(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Hello World (example publisher)

Description: This tutorial shows step by step how to create a publisher using rosserial.

Keywords: MBED, rosserial, serial

Tutorial Level: BEGINNER

Next Tutorial: Blink (example subscriber)

  Show EOL distros: 

Hello World: Creating a Publisher

The Code

We'll start our exploration into rosserial by creating a "hello world" program for our MBED. It is included as part of the examples for the MBED plataform of the rosserial repository.

Open the Hello World example placed on your previously downloaded rosserial/rosserial_mbed/examples directory, and open the HelloWorld.cpp file in your favorite text editor:

  •    1 /*
       2  * rosserial Publisher Example
       3  * Prints "hello world!"
       4  */
       5 
       6 #include"mbed.h"
       7 #include <ros.h>
       8 #include <std_msgs/String.h>
       9 
      10 ros::NodeHandle  nh;
      11 
      12 std_msgs::String str_msg;
      13 ros::Publisher chatter("chatter", &str_msg);
      14 
      15 char hello[13] = "hello world!";
      16 
      17 DigitalOut led = LED1;
      18 
      19 int main() {
      20     nh.initNode();
      21     nh.advertise(chatter);
      22 
      23     while (1) {
      24         led = !led;
      25         str_msg.data = hello;
      26         chatter.publish( &str_msg );
      27         nh.spinOnce();
      28         wait_ms(1000);
      29     }
      30 }
    

If you're using the official online compiler you can import this program using this link.

The Code Explained

Now, let's break the code down.

   6 #include"mbed.h"
   7 #include <ros.h>
   8 #include <std_msgs/String.h>
   9 

As a part of every ROS MBED program, you need to include the ros.h header file and header files for any messages that you will be using.

  10 ros::NodeHandle  nh;

Next, we need to instantiate the node handle, which allows our program to create publishers and subscribers. The node handle also takes care of serial port communications.

  12 std_msgs::String str_msg;
  13 ros::Publisher chatter("chatter", &str_msg);

We need to instantiate the publishers and subscribers that we will be using. Here we instantiate a Publisher with a topic name of "chatter". The second parameter to Publisher is a reference to the message instance to be used for publishing.

  20     nh.initNode();
  21     nh.advertise(chatter);

We need to initialize your ROS node handle, advertise any topics being published, and subscribe to any topics you wish to listen to.

  23     while (1) {
  24         led = !led;
  25         str_msg.data = hello;
  26         chatter.publish( &str_msg );
  27         nh.spinOnce();
  28         wait_ms(1000);
  29     }

Finally, inside the main function there's a loop, the node publishes "Hello World" and calls ros::spinOnce() where all of the ROS communication callbacks are handled, also there's a LED switching its state for every loop cycle.

Compiling and uploading the Code

As seen on the previous tutorial, you must compile the source code by using the makefile in order to generate the .bin file that will be uploaded later to your MBED board. This is no different from uploading any other mbed binary.

Running the Code

Now, launch the roscore in a new terminal window:

  • $ roscore

Next, run the rosserial client application that forwards your MBED messages to the rest of ROS. Make sure to use the correct serial port:

  • $ rosrun rosserial_python serial_node.py /dev/ttyACM0

Finally, watch the greetings come in from your MBED by launching a new terminal window and entering :

  • $ rostopic echo chatter

Further Reading

Please see rosserial/Overview for more information on publishers and subscribers. Also see limitations for information about more complex data types.

Wiki: rosserial_mbed/Tutorials/Hello World (last edited 2016-04-19 21:39:23 by GaryServin)